(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Getting Started with teer

Description: This tutorial guides you through the very first steps of using teer.

Tutorial Level: BEGINNER

Next Tutorial: Multiple Tasks

Why learn teer?

Teer, which stands for task-execution environment for robotics, is a Python library proposing the use of co-routines (called tasks) to implement executives. Teer is an alternative to executives based on state machines such as smach. Teer provides the following features:

  • Tasks are written as sequential code in standard Python.
  • Tasks can wait for a certain duration, for conditions to become true or for the termination of other tasks.
  • Tasks can create new tasks and kill other tasks.
  • Tasks can pause or resume other tasks.
  • Tasks are implemented as continuations (co-routines) using the Python yield keyword.

  • Conditions are evaluated as rarely as possible, avoiding regular polling of their expressions.
  • Waits use rospy.Time and rospy.Timer.

Compared to state-machines, teer allows to maintain sequential code for sequential actions, using multiple lightweight tasks to implement parallel flows of execution. Compared to multi-threading, the cooperative aspect of co-routines removes synchronisation hazards.

How to get more information

You can read the documentation on this wiki and the docstring. If you still have a question, you can ask it on answers.ros.org.

Creating your first task

Let us create our first task. Create a Python package as explained in the creating-package tutorial and put teer_ros, roslib and rospy as dependency. Call your package teer_tutorials and create a file named nodes/teer_getting_started.py in it. The first thing you have to do is to import the libraries:

   1 #!/usr/bin/env python
   2 import roslib; roslib.load_manifest('teer_tutorials')
   3 import rospy
   4 from teer_ros import *

A task in teer is a continuation, that is, a representation of the control state of a program. When you create a task, you have to give it a function that will be executed in the task's context. Before creating a task, you need to instantiate a Scheduler. The scheduler is responsible for managing tasks and running them. Let us create a scheduler and a function called hello_world(). For a function to be usable in a task, it must call yield at least one, to give the hand to the scheduler. If it does not, then there is no reason for it to be a task and not a normal function. To create a task, call the new_task function on the scheduler. This function returns the task identifier, which is the number you use to refer to the task when talking with scheduler:

   1 def hello_world():
   2     yield Pass()
   3     print('hello world!')
   4 
   5 rospy.init_node('teer_getting_started')
   6 sched = Scheduler()
   7 sched.new_task(hello_world())
   8 sched.run()

You should see that a task has been created, then hello world! printed, and then that the task has been terminated.

This task is not particularly interesting, so imagine that you want to wait 5 seconds between hello and world, you can change hello_world() to:

   1 def hello_world():
   2     print('hello')
   3     yield WaitDuration(5)
   4     print('world!')

You should see a wait of 5 seconds between hello and world. During this time, the task was suspended and the scheduler could run other tasks. We will see how to run multiple tasks in the next tutorial.

Wiki: executive_teer/Tutorials/Getting Started (last edited 2012-02-24 14:07:09 by StephaneMagnenat)